Class YoloObjectDetector

Class Documentation

class YoloObjectDetector

The core class for multiple object classification, detection and tracking.

Public Functions

explicit YoloObjectDetector()

Constructor.

~YoloObjectDetector()

Destructor. Free the reserved GPU memory.

void cameraCallback(const sensor_msgs::ImageConstPtr &image1, const sensor_msgs::ImageConstPtr &image2)

Callback for camera images published in ROS. In this function the ROS image ROS messages for left anf right view are stored in to OpenCV cv::Mat container and pad the images to be divisible by 4 to support stereo matching.

Parameters
  • image1 – Left image ROS message

  • image2 – Right image ROS message

cv::Mat getDepth(cv::Mat &leftFrame, cv::Mat &rightFrame)

This function returns the disparity image calculated using SGBM (Semi Global Block Matching) stereo matching algorithm.

Parameters
  • leftFrame – Rectified left camera view in grayscale. Image should be CV_8UC1 format. Width anf height of the image should be divisible by 4.

  • rightFrame – Rectified right camera view in grayscale. Image should be CV_8UC1 format. Width anf height of the image should be divisible by 4.

Returns

Disparity image in CV_8UC1 format. Disparity values are in the range of 0 to ‘disp_size’ (Defined in demo.launch under argument name ‘disparity_scope’, should either be 64 or 128).

void loadCameraCalibration(const sensor_msgs::CameraInfoConstPtr &left_info, const sensor_msgs::CameraInfoConstPtr &right_info)

In this function external and internal stereo camera parameters are read from ROS messages. ObstacleDetector class which is used to calculate obstacle points, road and slope is initialized.

Parameters
  • left_info – ROS message containing information on left camera and left images

  • right_info – ROS message containing information on right camera and right images

void DefineLUTs()

This function defines look up tables that stores 3D information (Z_depth, X_direction, Y_direction) for all the possible points and disparities for the quick access.

bool readParameters(ros::NodeHandle nh, ros::NodeHandle nh_p)

Reads and verifies the ROS parameters and parameters required for this code. (Parameters can be set in ‘demo.launch’ file)

Returns

true if successful.

Public Members

cv::Mat disparityFrame

Contains the current disparity image of type cv::Mat CV_8UC1. This is used in many functions when 3D information is required.

int globalframe
int Scale

This parameter is used to scale down the calibration parameters and image size and is a user input in the demo.launch file.

double stereo_baseline_

Baseline of the stereo rig.

double u0

Camera center in x-direction in the rectified image coordinates.

double v0

Camera center in y-direction in the rectified image coordinates.

double focal

Focal length of the rectified stereo rig.